[Documentation] [TitleIndex] [WordIndex

Only released in EOL distros:  

Package Summary

Dynamixel and 3mxl driver

Package Summary

Dynamixel and 3mxl driver

Documentation

Driver for Dynamixel servos and 3mxl motor board. This package provides a library and interactive test node, no ROS interface.

For the main API, see the documentation of the C3mxl class.

Initialization

Direct communication

You can either communicate using the standard Linux serial port API (/dev/ttyXXXX) or directly using the FTDI driver (if you have an FTDI USB to serial converter). The latter is generally faster and more reliable.

LxSerial

   1 #include <threemxl/C3mxl.h>
   2 
   3 // ...
   4 
   5 C3mxl *motor = new C3mxl();
   6 LxSerial *serial_port = new LxSerial();
   7 CDxlConfig *config = new CDxlConfig();
   8 
   9 serial_port->port_open("/dev/ttyUSB0", LxSerial::RS485_FTDI);
  10 serial_port->set_speed(LxSerial::S921600);
  11 motor->setSerialPort(serial_port);
  12 
  13 motor->setConfig(config->setID(109));
  14 motor->init(false);

LxFTDI

You can find the USB ID using lsusb.

   1 #include <threemxl/C3mxl.h>
   2 #include <threemxl/LxFTDI.h>
   3 
   4 // ...
   5 
   6 C3mxl *motor = new C3mxl();
   7 LxSerial *serial_port = new LxFTDI();
   8 CDxlConfig *config = new CDxlConfig();
   9 
  10 serial_port->port_open("i:0x0403:0x6001", LxSerial::RS485_FTDI);
  11 serial_port->set_speed_int(921600);
  12 motor->setSerialPort(serial_port);
  13 
  14 motor->setConfig(config->setID(109));
  15 motor->init(false);

shared_serial

To use multiple 3mxl boards on a single bus, use the shared_serial node and C3mxlROS class. A launch file would look like this:

<launch>
        <node name="threemxl_com" pkg="shared_serial" type="server" output="screen">
                <param name="port_name" value="/dev/ttyUSB1"/>
                <param name="port_type" value="RS485_FTDI"/>
                <param name="baud_rate" value="921600"/>
        </node>
        <node name="dxl_ros_example" pkg="threemxl" type="example" args="threemxl_com" output="screen"/>
</launch>

The motor can then be initialized using

   1 #include <threemxl/C3mxlROS.h>
   2 
   3 // ...
   4 
   5 C3mxlROS *motor = new C3mxlROS("/threemxl_com");
   6 CDxlConfig *config = new CDxlConfig();
   7 
   8 motor->setConfig(config->setID(109));
   9 motor->init(false);

Reading state

For efficiency reasons, reading state information is split in two sets of functions, get...() and present...(). get...() functions retrieve the state from the motor, while present...() functions return the information to the caller. An example:

   1 ros::Rate loop_rate(10);
   2 motor->setPos(0);
   3 do
   4 {
   5   loop_rate.sleep();
   6   motor->getPos();
   7 } while (ros::ok() && fabs(motor->presentPos()) > 0.01);

It is possible to retrieve more than one piece of state information at the same time, e.g. using getState().

Frequently Asked Questions


2023-10-28 13:07