Dynamixel_driver

This package handles dynamixel motors communication through dynamixel sdk.
It provides an interface to dynamixel_sdk.

Dynamixel Driver Node

The ROS Node is made to:
  • Send commands to dynamixel motors
  • Receive dynamixel motors data

Parameters - Dynamixel Driver

Dynamixel Driver’s Parameters
Name Description
dxl_hardware_control_loop_frequency
control loop frequency.
Default: ‘100.0’
dxl_hardware_write_frequency
Write frequency.
Default: ‘50.0’
dxl_hardware_read_data_frequency
Read frequency.
Default: ‘15.0’
dxl_hardware_read_status_frequency
Read dynamixels status frequency.
Default: ‘0.5’
dxl_hardware_check_connection_frequency
Check dynamixels connection frequency.
Default: ‘2.0’
dxl_motor_id_list
list of dynamixels ID
Default: ‘[2,3,6]’
dxl_motor_type_list
list of dynamixels type
Default: ‘[“xl430”,”xl430”,”xl320”]’

Services - Dynamixel Driver

Dynamixel Driver Package Services
Name Message Type Description
niryo_robot/dynamixel_driver/set_dxl_leds SetInt Control dynamixel LED
niryo_robot/dynamixel_driver/send_custom_dxl_value dynamixel_driver/SendCustomDxlValue Send a custom dynamixel command

Dependencies - Dynamixel Driver

Services & Messages files - Dynamixel Driver

SendCustomDxlValue (Service)

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

int8 motor_type # 3 (XL-320) or 2 (XL-430)
uint8 id
int32 value
int32 reg_address
int32 byte_number
---
int32 status
string message

DxlMotorHardwareStatus (Message)

niryo_robot_msgs/MotorHeader motor_identity

uint32 temperature
float64 voltage
uint32 error
string error_msg

DxlMotorCommand (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

DxlArrayMotorHardwareStatus (Message)

std_msgs/Header header
dynamixel_driver/DxlMotorHardwareStatus[] motors_hw_status