TTL Driver

This package handles motors which communicate via the protocol TTL.
This package is based on the DXL SDK. It provides an interface to dynamixel_sdk.

TTL Driver Node (For only the development and debugging propose)

The ROS Node is made to:
  • Initialize TTL Interface.
  • Get configuration of motors and add to TTL Interface.

TTL Interface Core

It is instantiated in Niryo Robot Hardware Interface package.

It has been conceived to:
  • Initialize the TTL Interface (Interface used by other packages) and physical bus with the configurations.
  • Add, remove and monitor devices.
  • Start getting data and sending data on the physical bus.
  • Start ROS stuffs like services, topics.

It belongs to the ROS namespace: /niryo_robot/ttl_driver/.

Parameters - TTL Driver

Note

These configuration parameters are chosen and tested many times to work correctly. Please make sure that you understand what you do before editing these files.

TTL Driver’s Parameters
Name Description
ttl_hardware_control_loop_frequency
Frequency of the bus control loop.
Default: ‘240.0’
ttl_hardware_write_frequency
Writes frequency on the bus.
Default: ‘120.0’
ttl_hardware_read_data_frequency
Reads frequency on the bus.
Default: ‘120.0’
ttl_hardware_read_status_frequency
Reads frequency for device status on the bus.
Default: ‘0.7’
ttl_hardware_read_end_effector_frequency
Read frequency for End Effector’s status.
Default: ‘13.0’
bus_params/Baudrate
Baudrates of TTL bus
Default: ‘1000000’
bus_params/uart_device_name
Name of UART port using
Default: ‘/dev/ttyAMA0’

Dependencies - TTL Driver

Services - TTL Driver

TTL Driver Package Services
Name Message Type Description
niryo_robot/ttl_driver/set_dxl_leds SetInt Controls dynamixel LED
niryo_robot/ttl_driver/send_custom_value SendCustomValue Writes data at a custom register address of a given TTL device
niryo_robot/ttl_driver/read_custom_value ReadCustomValue Reads data at a custom register address of a given TTL device
niryo_robot/ttl_driver/read_pid_value ReadPIDValue Reads the PID of dxl motors
niryo_robot/ttl_driver/write_pid_value WritePIDValue Writes the PID for dxl motors
niryo_robot/ttl_driver/read_velocity_profile ReadVelocityProfile Reads velocity Profile for steppers
niryo_robot/ttl_driver/write_velocity_profile WriteVelocityProfile Writes velocity Profile for steppers

Services & Messages files - TTL Driver

SendCustomValue (Service)

# Check XL-320 and XL-430 reference doc for
# the complete register table

uint8 id
int32 value
int32 reg_address
int32 byte_number
---
int32 status
string message

ReadCustomValue (Service)

# Check XL-320 and XL-430 reference doc for
# the complete register table

uint8 id
int32 reg_address
int32 byte_number
---
int32 value
int32 status
string message

ReadPIDValue (Service)

# Check XL-XXX motors reference doc for
# the complete register table

uint8 id
---
uint16 pos_p_gain
uint16 pos_i_gain
uint16 pos_d_gain

uint16 vel_p_gain
uint16 vel_i_gain

uint16 ff1_gain
uint16 ff2_gain

int32 status
string message

WritePIDValue (Service)

# Check XL-XXX motors reference doc for
# the complete register table

uint8 id
---
uint16 pos_p_gain
uint16 pos_i_gain
uint16 pos_d_gain

uint16 vel_p_gain
uint16 vel_i_gain

uint16 ff1_gain
uint16 ff2_gain

int32 status
string message

ReadVelocityProfile (Service)

# Check stepper ttl reference doc for
# the complete register table

uint8 id
---
float64 v_start

float64 a_1
float64 v_1

float64 a_max
float64 v_max
float64 d_max

float64 d_1

float64 v_stop

int32 status
string message

WriteVelocityProfile (Service)

# Check stepper ttl reference doc for
# the complete register table

uint8 id

float64 v_start

float64 a_1
float64 v_1

float64 a_max
float64 v_max
float64 d_max

float64 d_1

float64 v_stop
---
int32 status
string message

MotorHardwareStatus (Message)

niryo_robot_msgs/MotorHeader motor_identity

string firmware_version
uint32 temperature
float64 voltage
uint32 error
string error_msg

MotorCommand (Message)

uint8 cmd_type
uint8 CMD_TYPE_POSITION=1
uint8 CMD_TYPE_VELOCITY=2
uint8 CMD_TYPE_EFFORT=3
uint8 CMD_TYPE_TORQUE=4

uint8[] motors_id
uint32[] params

ArrayMotorHardwareStatus (Message)

std_msgs/Header header
ttl_driver/MotorHardwareStatus[] motors_hw_status